Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

navigator: fix acceptance radius for multicopter #17661

Merged
merged 2 commits into from
Jun 2, 2021

Conversation

julianoes
Copy link
Contributor

This fixes a regression introduced in #16646 which meant that the acceptance radius was no longer used at all for multicopter, and instead only the NAV_ACC_RAD param was used.

With this change we use the acceptance radius of the mission item again if it is actually set (and not NAN) which we did not do before, and we only do that for multicopter.

Found while working on mavlink/MAVSDK#1443.

@julianoes julianoes requested review from dagar and sfuhrer May 27, 2021 08:57

// We use the acceptance radius of the mission item if it has been set (not NAN)
// but only for multicopter.
if (_navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can't this logic live inside of get_acceptance_radius()? We could again pass _mission_item.acceptance_radius as an argument.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I actually found the way it was before quite confusing. So get_acceptance_radius() had this overload but the overload was only used from this location, right?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Right. If one anyway only wants to take the acceptance radius from the param then using get_default_acceptance_radius() would be cleaner though no? And always pass _mission_item.acceptance_radius as argument of get_acceptance_radius()?

@dagar
Copy link
Member

dagar commented May 28, 2021

3/4 SITL tests failed in "Fly VTOL mission". They all seem like they completed, but never disarmed.
https://github.com/PX4/PX4-Autopilot/pull/17661/checks?check_run_id=2683283777
https://logs.px4.io/plot_app?log=fc21c152-75ab-486b-aa4c-c7e316567998

Screen Shot 2021-05-27 at 9 44 55 PM

Restarting to get more data.

@julianoes
Copy link
Contributor Author

I'll see if I can reproduce.

LorenzMeier
LorenzMeier previously approved these changes May 28, 2021

// We use the acceptance radius of the mission item if it has been set (not NAN)
// but only for multicopter.
if (_navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Right. If one anyway only wants to take the acceptance radius from the param then using get_default_acceptance_radius() would be cleaner though no? And always pass _mission_item.acceptance_radius as argument of get_acceptance_radius()?

// We use the acceptance radius of the mission item if it has been set (not NAN)
// but only for multicopter.
if (_navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING
&& PX4_ISFINITE(_mission_item.acceptance_radius) && _mission_item.acceptance_radius > 0.0f) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is a comparison >0.0f safer than >FLT_EPSILON?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Right, let me change that.

@LorenzMeier
Copy link
Member

@julianoes SITL tests continue to fail - is this a release blocker? It is not a core safety issue as we default to the param in many other places, but some use cases might rely on setting the acceptance radius manually.

@julianoes
Copy link
Contributor Author

@LorenzMeier it makes sense to get it in before the release and I think the CI error is unrelated:

MAVLink: critical: Preflight Fail: vertical velocity estimate not stable (system_impl.cpp:254)

This fixes a regression introduced in
#16646
which meant that the acceptance radius was no longer used at all for
multicopter, and instead only the NAV_ACC_RAD param was used.

With this change we use the acceptance radius of the mission item again
if it is actually set (and not NAN) which we did not do before, and we
only do that for multicopter.
This seems to slip in e.g. as part of the VTOL_LAND command.
@LorenzMeier LorenzMeier merged commit 1b67187 into master Jun 2, 2021
@LorenzMeier LorenzMeier deleted the pr-acceptance-radius branch June 2, 2021 05:28
@Kim-zhi-jiang
Copy link

Only my suggestion
VTOL need 3 ACC RAD 1 FC point way , 2 MC , 3 VTOL back start RAD, we only one NAV_ACC_RAD.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants